Real-time Performance and Trajectory Jitter Troubleshooting
Arm movements have noticeable hitches and jitter in real-time setup
Problem: When running MoveIt Pro drivers container in real-time on x86/Intel or ARM/Nvidia Jetson platforms, arm motions show noticeable hitches and jitter that can be seen and felt during movement, even with real-time kernel and priority settings configured.
Solution: This issue typically manifests in two different ways that require different solutions:
For Large Jerky Motions (Real-time Performance Issues)
If you see large, irregular jerky motions, this indicates real-time performance problems. Try these Docker container CPU optimization settings in your docker-compose.yaml
:
services:
drivers:
# ... existing configuration ...
# Ensures the drivers container has RT priority
ulimits:
rtprio: 99
# CPU optimization options
cpuset-cpus: "0-3" # Pin to specific CPUs for isolation
cpu-shares: 2048 # Increase CPU priority (>1024)
For advanced real-time optimization, consider CPU isolation using boot parameters:
# Add to boot parameters
isolcpus=0,1 nohz_full=0,1 rcu_nocbs=0,1
Then pin the drivers container to those isolated CPUs:
services:
drivers:
cpuset-cpus: "0,1" # Use isolated CPUs
For Small Regular "Staccato" Jitter (Trajectory Configuration Issues)
If you see small, regular jitter where the arm appears to go to zero velocity at each trajectory step (creating a staccato effect), this is likely a trajectory configuration issue, not a real-time performance problem.
This can be caused by using both position and velocity command interfaces simultaneously. To fix this:
- Remove the velocity
command_interface
from yourros_controllers.yaml
file - Remove the velocity
command_interface
from your robot'sros2_control
xacro file - Ensure only the position command interface is used for joints
You can also try increasing the collision_check_rate
parameter in your MoveIt Servo YAML configuration to match your robot's duty cycle:
collision_check_rate: 100.0 # [Hz] Match your robot's expected duty cycle
If real-time optimization eliminates large jerky motions but small regular jitter persists, you've likely resolved the real-time issues and should focus on trajectory configuration instead.